(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Getting started with NXT leJOS, using nxt_lejos_proxy

Description: Getting started with NXT leJOS, using nxt_lejos_proxy

Keywords: NXT

Tutorial Level: BEGINNER

Installation

See nxt_lejos/Installation

Testing a Sensor

Before we start running a whole robot, let's take a first small step. Take your brick and attach an ultrasonic sensor to PORT 1.

Create a Scratch Package

Before starting this tutorial, take the time to create a scratch package to work in and manipulate the example code. See creating a ROS package to learn more about creating a package. In the nxt_lejos folder, create a package called learning_nxt_lejos, with a dependency on nxt_lejos_proxy:

  • roscd nxt_lejos
    roscreate-pkg learning_nxt_lejos nxt_lejos_proxy
    cd learning_nxt_lejos
    rm Makefile CMakeLists.txt

Configuration file

The nxt_lejos_proxy bindings need to know which sensors are connected to your brick, and which port they are connected to. This is described in a configuration file. For our example with only one sensor, let's create a configuration file called NXT.yaml that looks like this:

  • nxt_robot:
      - type: ultrasonic
        name: ultrasonic_sensor
        port: PORT_1
        desired_frequency: 20.0

This configuration tells nxt_lejos_proxy that we have on sensor which is an ultrasonic sensor. We give the sensor a name ultrasonic_sensor, and connect this sensor to PORT_1 on the brick. The desired frequency specifies how many times per second (Hz) we want to read the status of the ultrasonic sensor. Note that you can't set this frequency to some really big number, because the brick can't handle really high frequencies. 10 - 60Hz is typically a good value.

Launch file

Now all we need to do is create a ROS launch file that will start up nxt_lejos_ros. Let's create a launch file called proxy.launch:

  • <launch>
    <rosparam command="load" file="$(find learning_nxt_lejos)/NXT.yaml" />
    <param name="brick_name" value="NOISY"/>
    <param name="connection" value="bluetooth"/>
    <node pkg="nxt_lejos_proxy" 
            type="nxt_lejos_proxy" 
            args="org.lejos.ros.nodes.ROSProxy" 
            name="nxt_lejos_proxy" 
            output="screen">        
    </node>    
    </launch>

Running the ROS Responder

You must run the leJOS sample, ROSResponder, on your NXT. Upload the sample to the NXT and make it the default program. After you switch on the NXT brick, press enter to run the default program, and ROSResponder will run.

Running the test

Now we are ready to run the test. First, turn on your brick, and the run:

  • roslaunch proxy.launch

You should see some output like this:

  • started roslaunch server http://localhost:60631/
    
    SUMMARY
    ========
    
    PARAMETERS
     * /rosversion
     * /connection
     * /rosdistro
     * /nxt_robot
     * /brick_name
    
    NODES
      /
        nxt_lejos_proxy (nxt_lejos_proxy/nxt_lejos_proxy)
    
    auto-starting new master
    
    process[master]: started with pid [11282]
    ROS_MASTER_URI=http://localhost:11311
    
    setting /run_id to 8cb6fafe-d7da-11e1-b791-001676aada6c
    process[rosout-1]: started with pid [11295]
    started core service [/rosout]
    process[nxt_lejos_proxy-2]: started with pid [11298]
    Loading node class: org.lejos.ros.nodes.ROSProxy
    27-Jul-2012 12:02:27 org.ros.internal.node.client.Registrar <init>
    INFO: MasterXmlRpcEndpoint URI: http://localhost:11311
    27-Jul-2012 12:02:27 org.ros.internal.node.client.Registrar onPublisherAdded
    INFO: Registering publisher: Publisher<PublisherDefinition<PublisherIdentifier<NodeIdentifier</nxt_lejos_proxy, http://localhost:56303/>, TopicIdentifier</rosout>>, Topic<TopicIdentifier</rosout>, TopicDescription<rosgraph_msgs/Log, acffd30cd6b6de30f120938c17c593fb>>>>
    27-Jul-2012 12:02:27 org.ros.internal.node.client.Registrar callMaster
    INFO: Response<Success, Registered [/nxt_lejos_proxy] as publisher of [/rosout], [http://localhost:55158/]>
    27-Jul-2012 12:02:27 org.ros.internal.node.topic.DefaultPublisher$1 onMasterRegistrationSuccess
    INFO: Publisher registered: Publisher<PublisherDefinition<PublisherIdentifier<NodeIdentifier</nxt_lejos_proxy, http://localhost:56303/>, TopicIdentifier</rosout>>, Topic<TopicIdentifier</rosout>, TopicDescription<rosgraph_msgs/Log, acffd30cd6b6de30f120938c17c593fb>>>>
    Brick name is NOISY
    Connection is bluetooth
    * Connecting with a NXT brick
    BlueCove version 2.1.0 on bluez
    ROS node connected to NXT brick NOISY
    Type is ultrasonic
    Name is ultrasonic_sensor
    Port is PORT_1
    Desired frequency is 20.0
    27-Jul-2012 12:02:30 org.ros.internal.node.client.Registrar onPublisherAdded
    INFO: Registering publisher: Publisher<PublisherDefinition<PublisherIdentifier<NodeIdentifier</nxt_lejos_proxy, http://localhost:56303/>, TopicIdentifier</ultrasonic_sensor>>, Topic<TopicIdentifier</ultrasonic_sensor>, TopicDescription<sensor_msgs/Range, c005c34273dc426c67a020a87bc24148>>>>
    27-Jul-2012 12:02:30 org.ros.internal.node.client.Registrar callMaster
    INFO: Response<Success, Registered [/nxt_lejos_proxy] as publisher of [/ultrasonic_sensor], []>
    27-Jul-2012 12:02:30 org.ros.internal.node.topic.DefaultPublisher$1 onMasterRegistrationSuccess
    INFO: Publisher registered: Publisher<PublisherDefinition<PublisherIdentifier<NodeIdentifier</nxt_lejos_proxy, http://localhost:56303/>, TopicIdentifier</ultrasonic_sensor>>, Topic<TopicIdentifier</ultrasonic_sensor>, TopicDescription<sensor_msgs/Range, c005c34273dc426c67a020a87bc24148>>>>
    27-Jul-2012 12:02:30 org.ros.internal.node.client.Registrar onSubscriberAdded
    INFO: Registering subscriber: Subscriber<Topic<TopicIdentifier</play_tone>, TopicDescription<nxt_lejos_msgs/Tone, e1d9b86aeb1932bcd48bbf7f748a6c8d>>>
    27-Jul-2012 12:02:30 org.ros.internal.node.client.Registrar callMaster
    INFO: Response<Success, Subscribed to [/play_tone], []>
    27-Jul-2012 12:02:30 org.ros.internal.node.topic.DefaultSubscriber$1 onMasterRegistrationSuccess
    INFO: Subscriber registered: Subscriber<Topic<TopicIdentifier</play_tone>, TopicDescription<nxt_lejos_msgs/Tone, e1d9b86aeb1932bcd48bbf7f748a6c8d>>>
    27-Jul-2012 12:02:30 org.ros.internal.node.client.Registrar onPublisherAdded
    INFO: Registering publisher: Publisher<PublisherDefinition<PublisherIdentifier<NodeIdentifier</nxt_lejos_proxy, http://localhost:56303/>, TopicIdentifier</battery>>, Topic<TopicIdentifier</battery>, TopicDescription<nxt_lejos_msgs/Battery, cd1e97d74e6d797b46bc5a51e820e6ae>>>>
    27-Jul-2012 12:02:30 org.ros.internal.node.client.Registrar callMaster
    INFO: Response<Success, Registered [/nxt_lejos_proxy] as publisher of [/battery], []>
    27-Jul-2012 12:02:30 org.ros.internal.node.topic.DefaultPublisher$1 onMasterRegistrationSuccess
    INFO: Publisher registered: Publisher<PublisherDefinition<PublisherIdentifier<NodeIdentifier</nxt_lejos_proxy, http://localhost:56303/>, TopicIdentifier</battery>>, Topic<TopicIdentifier</battery>, TopicDescription<nxt_lejos_msgs/Battery, cd1e97d74e6d797b46bc5a51e820e6ae>>>>

Seeing the sensor values

Now, you can see that the sensor is visible in ROS. Type in a new terminal

  • rostopic list

You can see that ultrasonic_sensor is in the list!

To get the output of the touch sensor, run:

  • rostopic echo ultrasonic_sensor

Move the ultrasonic sensor around and point it at obstacles. See the range value change.

Wiki: nxt_lejos_proxy/Tutorials/Getting Started (last edited 2012-07-27 11:27:37 by LawrieGriffiths)